diff --git a/mavlink_lib/gemini/gemini.h b/mavlink_lib/gemini/gemini.h index 289076da6a4250f5436d00ebe66e1761a22aab68..af702ed5cb0c43f2ef1f0a0ef154a68b88605c98 100644 --- a/mavlink_lib/gemini/gemini.h +++ b/mavlink_lib/gemini/gemini.h @@ -11,7 +11,7 @@ #endif #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -186839194089598031 +#define MAVLINK_THIS_XML_HASH 5773125515893874178 #ifdef __cplusplus extern "C" { @@ -20,11 +20,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 9, 171, 162, 92, 76, 38, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_LENGTHS {0, 8, 1, 1, 1, 1, 5, 1, 1, 4, 4, 12, 8, 2, 4, 8, 1, 5, 5, 7, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 74, 64, 32, 44, 32, 32, 32, 32, 56, 21, 5, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 46, 28, 27, 53, 77, 9, 171, 162, 92, 76, 39, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 109, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 122, 141, 6, 245, 115, 43, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_CRCS {0, 136, 198, 165, 248, 184, 215, 160, 226, 113, 38, 71, 67, 218, 44, 81, 181, 110, 22, 65, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 50, 146, 57, 72, 87, 223, 245, 212, 140, 148, 6, 155, 87, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 109, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 242, 142, 108, 133, 234, 66, 122, 141, 6, 245, 115, 74, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} #endif #include "../protocol.h" @@ -180,6 +180,7 @@ typedef enum PinsList #include "./mavlink_msg_set_atomic_valve_timing_tc.h" #include "./mavlink_msg_set_valve_maximum_aperture_tc.h" #include "./mavlink_msg_conrig_state_tc.h" +#include "./mavlink_msg_set_ignition_time_tc.h" #include "./mavlink_msg_ack_tm.h" #include "./mavlink_msg_nack_tm.h" #include "./mavlink_msg_gps_tm.h" @@ -214,11 +215,11 @@ typedef enum PinsList #undef MAVLINK_THIS_XML_HASH -#define MAVLINK_THIS_XML_HASH -186839194089598031 +#define MAVLINK_THIS_XML_HASH 5773125515893874178 #if MAVLINK_THIS_XML_HASH == MAVLINK_PRIMARY_XML_HASH -# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_TARS_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TARS_TM", 207 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }} +# define MAVLINK_MESSAGE_INFO {{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING_TC, MAVLINK_MESSAGE_INFO_COMMAND_TC, MAVLINK_MESSAGE_INFO_SYSTEM_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SENSOR_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SERVO_TM_REQUEST_TC, MAVLINK_MESSAGE_INFO_SET_SERVO_ANGLE_TC, MAVLINK_MESSAGE_INFO_WIGGLE_SERVO_TC, MAVLINK_MESSAGE_INFO_RESET_SERVO_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_REFERENCE_TEMPERATURE_TC, MAVLINK_MESSAGE_INFO_SET_ORIENTATION_TC, MAVLINK_MESSAGE_INFO_SET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_RAW_EVENT_TC, MAVLINK_MESSAGE_INFO_SET_DEPLOYMENT_ALTITUDE_TC, MAVLINK_MESSAGE_INFO_SET_TARGET_COORDINATES_TC, MAVLINK_MESSAGE_INFO_SET_ALGORITHM_TC, MAVLINK_MESSAGE_INFO_SET_ATOMIC_VALVE_TIMING_TC, MAVLINK_MESSAGE_INFO_SET_VALVE_MAXIMUM_APERTURE_TC, MAVLINK_MESSAGE_INFO_CONRIG_STATE_TC, MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACK_TM, MAVLINK_MESSAGE_INFO_NACK_TM, MAVLINK_MESSAGE_INFO_GPS_TM, MAVLINK_MESSAGE_INFO_IMU_TM, MAVLINK_MESSAGE_INFO_PRESSURE_TM, MAVLINK_MESSAGE_INFO_ADC_TM, MAVLINK_MESSAGE_INFO_VOLTAGE_TM, MAVLINK_MESSAGE_INFO_CURRENT_TM, MAVLINK_MESSAGE_INFO_TEMP_TM, MAVLINK_MESSAGE_INFO_LOAD_TM, MAVLINK_MESSAGE_INFO_ATTITUDE_TM, MAVLINK_MESSAGE_INFO_SENSOR_STATE_TM, MAVLINK_MESSAGE_INFO_SERVO_TM, MAVLINK_MESSAGE_INFO_PIN_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_RECEIVER_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_TM, MAVLINK_MESSAGE_INFO_FSM_TM, MAVLINK_MESSAGE_INFO_LOGGER_TM, MAVLINK_MESSAGE_INFO_MAVLINK_STATS_TM, MAVLINK_MESSAGE_INFO_TASK_STATS_TM, MAVLINK_MESSAGE_INFO_ADA_TM, MAVLINK_MESSAGE_INFO_NAS_TM, MAVLINK_MESSAGE_INFO_TARS_TM, MAVLINK_MESSAGE_INFO_ROCKET_FLIGHT_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_FLIGHT_TM, MAVLINK_MESSAGE_INFO_ROCKET_STATS_TM, MAVLINK_MESSAGE_INFO_PAYLOAD_STATS_TM, MAVLINK_MESSAGE_INFO_GSE_TM, MAVLINK_MESSAGE_INFO_MOTOR_TM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +# define MAVLINK_MESSAGE_NAMES {{ "ACK_TM", 100 }, { "ADA_TM", 205 }, { "ADC_TM", 105 }, { "ATTITUDE_TM", 110 }, { "COMMAND_TC", 2 }, { "CONRIG_STATE_TC", 19 }, { "CURRENT_TM", 107 }, { "FSM_TM", 201 }, { "GPS_TM", 102 }, { "GSE_TM", 212 }, { "IMU_TM", 103 }, { "LOAD_TM", 109 }, { "LOGGER_TM", 202 }, { "MAVLINK_STATS_TM", 203 }, { "MOTOR_TM", 213 }, { "NACK_TM", 101 }, { "NAS_TM", 206 }, { "PAYLOAD_FLIGHT_TM", 209 }, { "PAYLOAD_STATS_TM", 211 }, { "PING_TC", 1 }, { "PIN_TM", 113 }, { "PRESSURE_TM", 104 }, { "RAW_EVENT_TC", 13 }, { "RECEIVER_TM", 150 }, { "RESET_SERVO_TC", 8 }, { "ROCKET_FLIGHT_TM", 208 }, { "ROCKET_STATS_TM", 210 }, { "SENSOR_STATE_TM", 111 }, { "SENSOR_TM_REQUEST_TC", 4 }, { "SERVO_TM", 112 }, { "SERVO_TM_REQUEST_TC", 5 }, { "SET_ALGORITHM_TC", 16 }, { "SET_ATOMIC_VALVE_TIMING_TC", 17 }, { "SET_COORDINATES_TC", 12 }, { "SET_DEPLOYMENT_ALTITUDE_TC", 14 }, { "SET_IGNITION_TIME_TC", 20 }, { "SET_ORIENTATION_TC", 11 }, { "SET_REFERENCE_ALTITUDE_TC", 9 }, { "SET_REFERENCE_TEMPERATURE_TC", 10 }, { "SET_SERVO_ANGLE_TC", 6 }, { "SET_TARGET_COORDINATES_TC", 15 }, { "SET_VALVE_MAXIMUM_APERTURE_TC", 18 }, { "SYSTEM_TM_REQUEST_TC", 3 }, { "SYS_TM", 200 }, { "TARS_TM", 207 }, { "TASK_STATS_TM", 204 }, { "TEMP_TM", 108 }, { "VOLTAGE_TM", 106 }, { "WIGGLE_SERVO_TC", 7 }} # if MAVLINK_COMMAND_24BIT # include "../mavlink_get_info.h" # endif diff --git a/mavlink_lib/gemini/mavlink.h b/mavlink_lib/gemini/mavlink.h index aac8dec9e53e3a1a91097377766663d3e9be5f06..01d41a64efea70d33aec6464319ec6772eed3b37 100644 --- a/mavlink_lib/gemini/mavlink.h +++ b/mavlink_lib/gemini/mavlink.h @@ -6,7 +6,7 @@ #ifndef MAVLINK_H #define MAVLINK_H -#define MAVLINK_PRIMARY_XML_HASH -186839194089598031 +#define MAVLINK_PRIMARY_XML_HASH 5773125515893874178 #ifndef MAVLINK_STX #define MAVLINK_STX 254 diff --git a/mavlink_lib/gemini/mavlink_msg_gse_tm.h b/mavlink_lib/gemini/mavlink_msg_gse_tm.h index 13987102f391bfafaa8b3ec215897cef816910e1..a9ebf4f261b7a91844cf937a968181ef15e686fe 100644 --- a/mavlink_lib/gemini/mavlink_msg_gse_tm.h +++ b/mavlink_lib/gemini/mavlink_msg_gse_tm.h @@ -15,18 +15,19 @@ typedef struct __mavlink_gse_tm_t { uint8_t arming_state; /*< 1 If the rocket is armed*/ uint8_t filling_valve_state; /*< 1 If the filling valve is open*/ uint8_t venting_valve_state; /*< 1 If the venting valve is open*/ - uint8_t release_vlave_state; /*< 1 If the release valve is open*/ + uint8_t release_valve_state; /*< 1 If the release valve is open*/ + uint8_t main_valve_state; /*< 1 If the main valve is open */ uint8_t ignition_state; /*< 1 If the RIG is in ignition process*/ uint8_t tars_state; /*< 1 If the TARS algorithm is running*/ } mavlink_gse_tm_t; -#define MAVLINK_MSG_ID_GSE_TM_LEN 38 -#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 38 -#define MAVLINK_MSG_ID_212_LEN 38 -#define MAVLINK_MSG_ID_212_MIN_LEN 38 +#define MAVLINK_MSG_ID_GSE_TM_LEN 39 +#define MAVLINK_MSG_ID_GSE_TM_MIN_LEN 39 +#define MAVLINK_MSG_ID_212_LEN 39 +#define MAVLINK_MSG_ID_212_MIN_LEN 39 -#define MAVLINK_MSG_ID_GSE_TM_CRC 43 -#define MAVLINK_MSG_ID_212_CRC 43 +#define MAVLINK_MSG_ID_GSE_TM_CRC 74 +#define MAVLINK_MSG_ID_212_CRC 74 @@ -34,7 +35,7 @@ typedef struct __mavlink_gse_tm_t { #define MAVLINK_MESSAGE_INFO_GSE_TM { \ 212, \ "GSE_TM", \ - 13, \ + 14, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \ { "loadcell_tank", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_tank) }, \ { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \ @@ -43,9 +44,10 @@ typedef struct __mavlink_gse_tm_t { { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \ { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \ { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \ - { "release_vlave_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_vlave_state) }, \ - { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, ignition_state) }, \ - { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, tars_state) }, \ + { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \ + { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \ + { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \ + { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \ { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \ { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \ } \ @@ -53,7 +55,7 @@ typedef struct __mavlink_gse_tm_t { #else #define MAVLINK_MESSAGE_INFO_GSE_TM { \ "GSE_TM", \ - 13, \ + 14, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gse_tm_t, timestamp) }, \ { "loadcell_tank", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gse_tm_t, loadcell_tank) }, \ { "loadcell_vessel", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gse_tm_t, loadcell_vessel) }, \ @@ -62,9 +64,10 @@ typedef struct __mavlink_gse_tm_t { { "arming_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gse_tm_t, arming_state) }, \ { "filling_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gse_tm_t, filling_valve_state) }, \ { "venting_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gse_tm_t, venting_valve_state) }, \ - { "release_vlave_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_vlave_state) }, \ - { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, ignition_state) }, \ - { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, tars_state) }, \ + { "release_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_gse_tm_t, release_valve_state) }, \ + { "main_valve_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gse_tm_t, main_valve_state) }, \ + { "ignition_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gse_tm_t, ignition_state) }, \ + { "tars_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gse_tm_t, tars_state) }, \ { "battery_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gse_tm_t, battery_voltage) }, \ { "current_consumption", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gse_tm_t, current_consumption) }, \ } \ @@ -85,7 +88,8 @@ typedef struct __mavlink_gse_tm_t { * @param arming_state 1 If the rocket is armed * @param filling_valve_state 1 If the filling valve is open * @param venting_valve_state 1 If the venting valve is open - * @param release_vlave_state 1 If the release valve is open + * @param release_valve_state 1 If the release valve is open + * @param main_valve_state 1 If the main valve is open * @param ignition_state 1 If the RIG is in ignition process * @param tars_state 1 If the TARS algorithm is running * @param battery_voltage Battery voltage @@ -93,7 +97,7 @@ typedef struct __mavlink_gse_tm_t { * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_vlave_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) + uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GSE_TM_LEN]; @@ -107,9 +111,10 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon _mav_put_uint8_t(buf, 32, arming_state); _mav_put_uint8_t(buf, 33, filling_valve_state); _mav_put_uint8_t(buf, 34, venting_valve_state); - _mav_put_uint8_t(buf, 35, release_vlave_state); - _mav_put_uint8_t(buf, 36, ignition_state); - _mav_put_uint8_t(buf, 37, tars_state); + _mav_put_uint8_t(buf, 35, release_valve_state); + _mav_put_uint8_t(buf, 36, main_valve_state); + _mav_put_uint8_t(buf, 37, ignition_state); + _mav_put_uint8_t(buf, 38, tars_state); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN); #else @@ -124,7 +129,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon packet.arming_state = arming_state; packet.filling_valve_state = filling_valve_state; packet.venting_valve_state = venting_valve_state; - packet.release_vlave_state = release_vlave_state; + packet.release_valve_state = release_valve_state; + packet.main_valve_state = main_valve_state; packet.ignition_state = ignition_state; packet.tars_state = tars_state; @@ -149,7 +155,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon * @param arming_state 1 If the rocket is armed * @param filling_valve_state 1 If the filling valve is open * @param venting_valve_state 1 If the venting valve is open - * @param release_vlave_state 1 If the release valve is open + * @param release_valve_state 1 If the release valve is open + * @param main_valve_state 1 If the main valve is open * @param ignition_state 1 If the RIG is in ignition process * @param tars_state 1 If the TARS algorithm is running * @param battery_voltage Battery voltage @@ -158,7 +165,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack(uint8_t system_id, uint8_t compon */ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t timestamp,float loadcell_tank,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_vlave_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption) + uint64_t timestamp,float loadcell_tank,float loadcell_vessel,float filling_pressure,float vessel_pressure,uint8_t arming_state,uint8_t filling_valve_state,uint8_t venting_valve_state,uint8_t release_valve_state,uint8_t main_valve_state,uint8_t ignition_state,uint8_t tars_state,float battery_voltage,float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GSE_TM_LEN]; @@ -172,9 +179,10 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c _mav_put_uint8_t(buf, 32, arming_state); _mav_put_uint8_t(buf, 33, filling_valve_state); _mav_put_uint8_t(buf, 34, venting_valve_state); - _mav_put_uint8_t(buf, 35, release_vlave_state); - _mav_put_uint8_t(buf, 36, ignition_state); - _mav_put_uint8_t(buf, 37, tars_state); + _mav_put_uint8_t(buf, 35, release_valve_state); + _mav_put_uint8_t(buf, 36, main_valve_state); + _mav_put_uint8_t(buf, 37, ignition_state); + _mav_put_uint8_t(buf, 38, tars_state); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GSE_TM_LEN); #else @@ -189,7 +197,8 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c packet.arming_state = arming_state; packet.filling_valve_state = filling_valve_state; packet.venting_valve_state = venting_valve_state; - packet.release_vlave_state = release_vlave_state; + packet.release_valve_state = release_valve_state; + packet.main_valve_state = main_valve_state; packet.ignition_state = ignition_state; packet.tars_state = tars_state; @@ -210,7 +219,7 @@ static inline uint16_t mavlink_msg_gse_tm_pack_chan(uint8_t system_id, uint8_t c */ static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm) { - return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_vlave_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); + return mavlink_msg_gse_tm_pack(system_id, component_id, msg, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); } /** @@ -224,7 +233,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode(uint8_t system_id, uint8_t comp */ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gse_tm_t* gse_tm) { - return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_vlave_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); + return mavlink_msg_gse_tm_pack_chan(system_id, component_id, chan, msg, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); } /** @@ -239,7 +248,8 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t * @param arming_state 1 If the rocket is armed * @param filling_valve_state 1 If the filling valve is open * @param venting_valve_state 1 If the venting valve is open - * @param release_vlave_state 1 If the release valve is open + * @param release_valve_state 1 If the release valve is open + * @param main_valve_state 1 If the main valve is open * @param ignition_state 1 If the RIG is in ignition process * @param tars_state 1 If the TARS algorithm is running * @param battery_voltage Battery voltage @@ -247,7 +257,7 @@ static inline uint16_t mavlink_msg_gse_tm_encode_chan(uint8_t system_id, uint8_t */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_vlave_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) +static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GSE_TM_LEN]; @@ -261,9 +271,10 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time _mav_put_uint8_t(buf, 32, arming_state); _mav_put_uint8_t(buf, 33, filling_valve_state); _mav_put_uint8_t(buf, 34, venting_valve_state); - _mav_put_uint8_t(buf, 35, release_vlave_state); - _mav_put_uint8_t(buf, 36, ignition_state); - _mav_put_uint8_t(buf, 37, tars_state); + _mav_put_uint8_t(buf, 35, release_valve_state); + _mav_put_uint8_t(buf, 36, main_valve_state); + _mav_put_uint8_t(buf, 37, ignition_state); + _mav_put_uint8_t(buf, 38, tars_state); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC); #else @@ -278,7 +289,8 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time packet.arming_state = arming_state; packet.filling_valve_state = filling_valve_state; packet.venting_valve_state = venting_valve_state; - packet.release_vlave_state = release_vlave_state; + packet.release_valve_state = release_valve_state; + packet.main_valve_state = main_valve_state; packet.ignition_state = ignition_state; packet.tars_state = tars_state; @@ -294,7 +306,7 @@ static inline void mavlink_msg_gse_tm_send(mavlink_channel_t chan, uint64_t time static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const mavlink_gse_tm_t* gse_tm) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_vlave_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); + mavlink_msg_gse_tm_send(chan, gse_tm->timestamp, gse_tm->loadcell_tank, gse_tm->loadcell_vessel, gse_tm->filling_pressure, gse_tm->vessel_pressure, gse_tm->arming_state, gse_tm->filling_valve_state, gse_tm->venting_valve_state, gse_tm->release_valve_state, gse_tm->main_valve_state, gse_tm->ignition_state, gse_tm->tars_state, gse_tm->battery_voltage, gse_tm->current_consumption); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, (const char *)gse_tm, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC); #endif @@ -308,7 +320,7 @@ static inline void mavlink_msg_gse_tm_send_struct(mavlink_channel_t chan, const is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_vlave_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) +static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float loadcell_tank, float loadcell_vessel, float filling_pressure, float vessel_pressure, uint8_t arming_state, uint8_t filling_valve_state, uint8_t venting_valve_state, uint8_t release_valve_state, uint8_t main_valve_state, uint8_t ignition_state, uint8_t tars_state, float battery_voltage, float current_consumption) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -322,9 +334,10 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin _mav_put_uint8_t(buf, 32, arming_state); _mav_put_uint8_t(buf, 33, filling_valve_state); _mav_put_uint8_t(buf, 34, venting_valve_state); - _mav_put_uint8_t(buf, 35, release_vlave_state); - _mav_put_uint8_t(buf, 36, ignition_state); - _mav_put_uint8_t(buf, 37, tars_state); + _mav_put_uint8_t(buf, 35, release_valve_state); + _mav_put_uint8_t(buf, 36, main_valve_state); + _mav_put_uint8_t(buf, 37, ignition_state); + _mav_put_uint8_t(buf, 38, tars_state); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GSE_TM, buf, MAVLINK_MSG_ID_GSE_TM_MIN_LEN, MAVLINK_MSG_ID_GSE_TM_LEN, MAVLINK_MSG_ID_GSE_TM_CRC); #else @@ -339,7 +352,8 @@ static inline void mavlink_msg_gse_tm_send_buf(mavlink_message_t *msgbuf, mavlin packet->arming_state = arming_state; packet->filling_valve_state = filling_valve_state; packet->venting_valve_state = venting_valve_state; - packet->release_vlave_state = release_vlave_state; + packet->release_valve_state = release_valve_state; + packet->main_valve_state = main_valve_state; packet->ignition_state = ignition_state; packet->tars_state = tars_state; @@ -434,15 +448,25 @@ static inline uint8_t mavlink_msg_gse_tm_get_venting_valve_state(const mavlink_m } /** - * @brief Get field release_vlave_state from gse_tm message + * @brief Get field release_valve_state from gse_tm message * * @return 1 If the release valve is open */ -static inline uint8_t mavlink_msg_gse_tm_get_release_vlave_state(const mavlink_message_t* msg) +static inline uint8_t mavlink_msg_gse_tm_get_release_valve_state(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 35); } +/** + * @brief Get field main_valve_state from gse_tm message + * + * @return 1 If the main valve is open + */ +static inline uint8_t mavlink_msg_gse_tm_get_main_valve_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + /** * @brief Get field ignition_state from gse_tm message * @@ -450,7 +474,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_release_vlave_state(const mavlink_m */ static inline uint8_t mavlink_msg_gse_tm_get_ignition_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 36); + return _MAV_RETURN_uint8_t(msg, 37); } /** @@ -460,7 +484,7 @@ static inline uint8_t mavlink_msg_gse_tm_get_ignition_state(const mavlink_messag */ static inline uint8_t mavlink_msg_gse_tm_get_tars_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 37); + return _MAV_RETURN_uint8_t(msg, 38); } /** @@ -502,7 +526,8 @@ static inline void mavlink_msg_gse_tm_decode(const mavlink_message_t* msg, mavli gse_tm->arming_state = mavlink_msg_gse_tm_get_arming_state(msg); gse_tm->filling_valve_state = mavlink_msg_gse_tm_get_filling_valve_state(msg); gse_tm->venting_valve_state = mavlink_msg_gse_tm_get_venting_valve_state(msg); - gse_tm->release_vlave_state = mavlink_msg_gse_tm_get_release_vlave_state(msg); + gse_tm->release_valve_state = mavlink_msg_gse_tm_get_release_valve_state(msg); + gse_tm->main_valve_state = mavlink_msg_gse_tm_get_main_valve_state(msg); gse_tm->ignition_state = mavlink_msg_gse_tm_get_ignition_state(msg); gse_tm->tars_state = mavlink_msg_gse_tm_get_tars_state(msg); #else diff --git a/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h b/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h index c668f830d94289c491a99441f44a0354bb6e54e5..767be290e5f5524ce02c1663f7eaedcd12a5a34f 100644 --- a/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h +++ b/mavlink_lib/gemini/mavlink_msg_set_atomic_valve_timing_tc.h @@ -5,7 +5,7 @@ typedef struct __mavlink_set_atomic_valve_timing_tc_t { - uint32_t maximum_timing; /*< Maximum timing in [sec]*/ + uint32_t maximum_timing; /*< [ms] Maximum timing in [ms]*/ uint8_t servo_id; /*< A member of the ServosList enum*/ } mavlink_set_atomic_valve_timing_tc_t; @@ -45,7 +45,7 @@ typedef struct __mavlink_set_atomic_valve_timing_tc_t { * @param msg The MAVLink message to compress the data into * * @param servo_id A member of the ServosList enum - * @param maximum_timing Maximum timing in [sec] + * @param maximum_timing [ms] Maximum timing in [ms] * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack(uint8_t syste * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param servo_id A member of the ServosList enum - * @param maximum_timing Maximum timing in [sec] + * @param maximum_timing [ms] Maximum timing in [ms] * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_set_atomic_valve_timing_tc_encode_chan(uint8_ * @param chan MAVLink channel to send the message * * @param servo_id A member of the ServosList enum - * @param maximum_timing Maximum timing in [sec] + * @param maximum_timing [ms] Maximum timing in [ms] */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -212,7 +212,7 @@ static inline uint8_t mavlink_msg_set_atomic_valve_timing_tc_get_servo_id(const /** * @brief Get field maximum_timing from set_atomic_valve_timing_tc message * - * @return Maximum timing in [sec] + * @return [ms] Maximum timing in [ms] */ static inline uint32_t mavlink_msg_set_atomic_valve_timing_tc_get_maximum_timing(const mavlink_message_t* msg) { diff --git a/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h b/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h new file mode 100644 index 0000000000000000000000000000000000000000..8ca91d61d9f9331adcf84943b20765cc5b65bc74 --- /dev/null +++ b/mavlink_lib/gemini/mavlink_msg_set_ignition_time_tc.h @@ -0,0 +1,213 @@ +#pragma once +// MESSAGE SET_IGNITION_TIME_TC PACKING + +#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC 20 + + +typedef struct __mavlink_set_ignition_time_tc_t { + uint32_t timing; /*< [ms] Timing in [ms]*/ +} mavlink_set_ignition_time_tc_t; + +#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN 4 +#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN 4 +#define MAVLINK_MSG_ID_20_LEN 4 +#define MAVLINK_MSG_ID_20_MIN_LEN 4 + +#define MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC 79 +#define MAVLINK_MSG_ID_20_CRC 79 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \ + 20, \ + "SET_IGNITION_TIME_TC", \ + 1, \ + { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_SET_IGNITION_TIME_TC { \ + "SET_IGNITION_TIME_TC", \ + 1, \ + { { "timing", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_ignition_time_tc_t, timing) }, \ + } \ +} +#endif + +/** + * @brief Pack a set_ignition_time_tc message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timing [ms] Timing in [ms] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_ignition_time_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t timing) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN]; + _mav_put_uint32_t(buf, 0, timing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN); +#else + mavlink_set_ignition_time_tc_t packet; + packet.timing = timing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +} + +/** + * @brief Pack a set_ignition_time_tc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timing [ms] Timing in [ms] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_ignition_time_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t timing) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN]; + _mav_put_uint32_t(buf, 0, timing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN); +#else + mavlink_set_ignition_time_tc_t packet; + packet.timing = timing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_IGNITION_TIME_TC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +} + +/** + * @brief Encode a set_ignition_time_tc struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_ignition_time_tc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_ignition_time_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc) +{ + return mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, msg, set_ignition_time_tc->timing); +} + +/** + * @brief Encode a set_ignition_time_tc struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_ignition_time_tc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_ignition_time_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc) +{ + return mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, chan, msg, set_ignition_time_tc->timing); +} + +/** + * @brief Send a set_ignition_time_tc message + * @param chan MAVLink channel to send the message + * + * @param timing [ms] Timing in [ms] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_ignition_time_tc_send(mavlink_channel_t chan, uint32_t timing) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN]; + _mav_put_uint32_t(buf, 0, timing); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +#else + mavlink_set_ignition_time_tc_t packet; + packet.timing = timing; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)&packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +#endif +} + +/** + * @brief Send a set_ignition_time_tc message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_set_ignition_time_tc_send_struct(mavlink_channel_t chan, const mavlink_set_ignition_time_tc_t* set_ignition_time_tc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_set_ignition_time_tc_send(chan, set_ignition_time_tc->timing); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)set_ignition_time_tc, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +#endif +} + +#if MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This variant of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_ignition_time_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timing) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, timing); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, buf, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +#else + mavlink_set_ignition_time_tc_t *packet = (mavlink_set_ignition_time_tc_t *)msgbuf; + packet->timing = timing; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC, (const char *)packet, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_CRC); +#endif +} +#endif + +#endif + +// MESSAGE SET_IGNITION_TIME_TC UNPACKING + + +/** + * @brief Get field timing from set_ignition_time_tc message + * + * @return [ms] Timing in [ms] + */ +static inline uint32_t mavlink_msg_set_ignition_time_tc_get_timing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a set_ignition_time_tc message into a struct + * + * @param msg The message to decode + * @param set_ignition_time_tc C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_ignition_time_tc_decode(const mavlink_message_t* msg, mavlink_set_ignition_time_tc_t* set_ignition_time_tc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + set_ignition_time_tc->timing = mavlink_msg_set_ignition_time_tc_get_timing(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN? msg->len : MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN; + memset(set_ignition_time_tc, 0, MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_LEN); + memcpy(set_ignition_time_tc, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/mavlink_lib/gemini/testsuite.h b/mavlink_lib/gemini/testsuite.h index e281f97153e3549b8798fd67ee1238574dfa6ce3..3a74cccc6004c94b7e0eab9c3fc0c4c788170196 100644 --- a/mavlink_lib/gemini/testsuite.h +++ b/mavlink_lib/gemini/testsuite.h @@ -1160,6 +1160,65 @@ static void mavlink_test_conrig_state_tc(uint8_t system_id, uint8_t component_id #endif } +static void mavlink_test_set_ignition_time_tc(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_SET_IGNITION_TIME_TC >= 256) { + return; + } +#endif + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_set_ignition_time_tc_t packet_in = { + 963497464 + }; + mavlink_set_ignition_time_tc_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.timing = packet_in.timing; + + +#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 + if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + // cope with extensions + memset(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_IGNITION_TIME_TC_MIN_LEN); + } +#endif + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_ignition_time_tc_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_ignition_time_tc_pack(system_id, component_id, &msg , packet1.timing ); + mavlink_msg_set_ignition_time_tc_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_ignition_time_tc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timing ); + mavlink_msg_set_ignition_time_tc_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_set_ignition_time_tc_decode(last_msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_ignition_time_tc_send(MAVLINK_COMM_1 , packet1.timing ); + mavlink_msg_set_ignition_time_tc_decode(last_msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + +#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO + MAVLINK_ASSERT(mavlink_get_message_info_by_name("SET_IGNITION_TIME_TC") != NULL); + MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_SET_IGNITION_TIME_TC) != NULL); +#endif +} + static void mavlink_test_ack_tm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) { #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 @@ -3015,7 +3074,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_gse_tm_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235,46,113,180 + 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,101,168,235,46,113,180,247 }; mavlink_gse_tm_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); @@ -3029,7 +3088,8 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink packet1.arming_state = packet_in.arming_state; packet1.filling_valve_state = packet_in.filling_valve_state; packet1.venting_valve_state = packet_in.venting_valve_state; - packet1.release_vlave_state = packet_in.release_vlave_state; + packet1.release_valve_state = packet_in.release_valve_state; + packet1.main_valve_state = packet_in.main_valve_state; packet1.ignition_state = packet_in.ignition_state; packet1.tars_state = packet_in.tars_state; @@ -3046,12 +3106,12 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_vlave_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); + mavlink_msg_gse_tm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_gse_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_vlave_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); + mavlink_msg_gse_tm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_gse_tm_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3064,7 +3124,7 @@ static void mavlink_test_gse_tm(uint8_t system_id, uint8_t component_id, mavlink MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_vlave_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); + mavlink_msg_gse_tm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.loadcell_tank , packet1.loadcell_vessel , packet1.filling_pressure , packet1.vessel_pressure , packet1.arming_state , packet1.filling_valve_state , packet1.venting_valve_state , packet1.release_valve_state , packet1.main_valve_state , packet1.ignition_state , packet1.tars_state , packet1.battery_voltage , packet1.current_consumption ); mavlink_msg_gse_tm_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3160,6 +3220,7 @@ static void mavlink_test_gemini(uint8_t system_id, uint8_t component_id, mavlink mavlink_test_set_atomic_valve_timing_tc(system_id, component_id, last_msg); mavlink_test_set_valve_maximum_aperture_tc(system_id, component_id, last_msg); mavlink_test_conrig_state_tc(system_id, component_id, last_msg); + mavlink_test_set_ignition_time_tc(system_id, component_id, last_msg); mavlink_test_ack_tm(system_id, component_id, last_msg); mavlink_test_nack_tm(system_id, component_id, last_msg); mavlink_test_gps_tm(system_id, component_id, last_msg); diff --git a/mavlink_lib/gemini/version.h b/mavlink_lib/gemini/version.h index 1fd61d311c9a9c71584a8814819875e22c3f5f02..60862b8d4c36fb6ce895b431c43cc05b5c3c6fb8 100644 --- a/mavlink_lib/gemini/version.h +++ b/mavlink_lib/gemini/version.h @@ -7,7 +7,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sat Apr 15 2023" +#define MAVLINK_BUILD_DATE "Fri Apr 21 2023" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 171 diff --git a/message_definitions/gemini.xml b/message_definitions/gemini.xml index 98513a6f6ff4062c41ad1ee59af089de06744fbf..8f5f27ee59d0e1daec1adea313720245ec0914d8 100644 --- a/message_definitions/gemini.xml +++ b/message_definitions/gemini.xml @@ -284,7 +284,7 @@ <message id="17" name="SET_ATOMIC_VALVE_TIMING_TC"> <description>Sets the maximum time that the valves can be open atomically</description> <field name="servo_id" type="uint8_t">A member of the ServosList enum</field> - <field name="maximum_timing" type="uint32_t">Maximum timing in [ms]</field> + <field name="maximum_timing" type="uint32_t" units="ms">Maximum timing in [ms]</field> </message> <message id="18" name="SET_VALVE_MAXIMUM_APERTURE_TC"> <description>Sets the maximum aperture of the specified valve. Set as value from 0 to 1</description> @@ -301,6 +301,10 @@ <field name="start_tars_btn" type="uint8_t">Startup TARS pressed</field> <field name="arm_switch" type="uint8_t">Arming switch state</field> </message> + <message id="20" name="SET_IGNITION_TIME_TC"> + <description>Sets the time in ms that the igniter stays on before the oxidant valve is opened</description> + <field name="timing" type="uint32_t" units="ms">Timing in [ms]</field> + </message> <!-- FROM ROCKET TO GROUND: GENERIC --> <message id="100" name="ACK_TM"> @@ -676,7 +680,8 @@ <field name="arming_state" type="uint8_t">1 If the rocket is armed</field> <field name="filling_valve_state" type="uint8_t">1 If the filling valve is open</field> <field name="venting_valve_state" type="uint8_t">1 If the venting valve is open</field> - <field name="release_vlave_state" type="uint8_t">1 If the release valve is open</field> + <field name="release_valve_state" type="uint8_t">1 If the release valve is open</field> + <field name="main_valve_state" type="uint8_t"> 1 If the main valve is open </field> <field name="ignition_state" type="uint8_t">1 If the RIG is in ignition process</field> <field name="tars_state" type="uint8_t">1 If the TARS algorithm is running</field> <field name="battery_voltage" type="float">Battery voltage</field>