diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 0575757a92..ce74664672 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1856,8 +1856,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) gcs[chan-MAVLINK_COMM_0].send_autopilot_version(); break; - case MAVLINK_MSG_ID_LED_CONTROL: - // send message to Notify + case MAVLINK_MSG_ID_LED_CONTROL_PATTERN: + case MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM: + case MAVLINK_MSG_ID_LED_CONTROL_MACRO: + // send message to AP_Notify AP_Notify::handle_led_control(msg); break; diff --git a/libraries/AP_Notify/OreoLED_PX4.cpp b/libraries/AP_Notify/OreoLED_PX4.cpp index 3b15f7657e..9386493c9c 100644 --- a/libraries/AP_Notify/OreoLED_PX4.cpp +++ b/libraries/AP_Notify/OreoLED_PX4.cpp @@ -45,11 +45,14 @@ OreoLED_PX4::OreoLED_PX4() : NotifyDevice(), _oreoled_fd(-1), _send_required(false), _state_desired_semaphore(false), - _pattern_override(0) + _mavlink_override(false) { // initialise desired and sent state memset(_state_desired,0,sizeof(_state_desired)); memset(_state_sent,0,sizeof(_state_sent)); + + memset(_desired_pattern, 0, sizeof(_desired_pattern)); + memset(_desired_param_update, 0, sizeof(_desired_param_update)); } // init - initialised the device @@ -91,14 +94,7 @@ void OreoLED_PX4::update() if (AP_Notify::flags.firmware_update) { // Force a syncronisation before setting the free-running colour cycle macro send_sync(); - set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_COLOUR_CYCLE); - return; - } - - // return immediately if custom pattern has been sent - if (OreoLED_PX4::_pattern_override != 0) { - // reset stage so patterns will be resent once override clears - last_stage = 0; + set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_FWUPDATE); return; } @@ -109,6 +105,13 @@ void OreoLED_PX4::update() } counter = 0; + // return immediately if custom pattern has been sent + if (_mavlink_override) { + // reset stage so patterns will be resent once override clears + last_stage = 0; + return; + } + // move forward one step step++; if (step >= 10) { @@ -207,7 +210,7 @@ void OreoLED_PX4::update() if (AP_Notify::flags.autopilot_mode) { // autopilot flight modes start breathing macro set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_AUTOMOBILE); - set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_BREATH); + set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_BREATHE); } else { // manual flight modes stop breathing -- solid color set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_AUTOMOBILE); @@ -220,6 +223,76 @@ void OreoLED_PX4::update() } } +// set_pattern - set a pattern with all parameters +void OreoLED_PX4::set_pattern(oreoled_patternset_t *pattern_args) +{ + // return immediately if no healty leds + if (!_overall_health) { + return; + } + + // get semaphore + _state_desired_semaphore = true; + + // check for all instances + if (pattern_args->instance == OREOLED_INSTANCE_ALL) { + // store desired pattern for all LEDs + for (uint8_t i = 0; i < OREOLED_NUM_LEDS; i++) { + if (_state_desired[i].mode != OREOLED_MODE_PATTERN) { + _state_desired[i].mode = OREOLED_MODE_PATTERN; + memcpy(&_desired_pattern[i], pattern_args, sizeof(_desired_pattern[0])); + _desired_pattern[i].instance = i; + } + } + _send_required = true; + } else if (pattern_args->instance < OREOLED_NUM_LEDS) { + // store desired pattern for one LED + if (_state_desired[pattern_args->instance].mode != OREOLED_MODE_PATTERN) { + _state_desired[pattern_args->instance].mode = OREOLED_MODE_PATTERN; + memcpy(&_desired_pattern[pattern_args->instance], pattern_args, sizeof(_desired_pattern[0])); + } + _send_required = true; + } + + // release semaphore + _state_desired_semaphore = false; +} + +// set_pattern_param - set an individual pattern parameter +void OreoLED_PX4::set_pattern_param(oreoled_paramupdate_t *paramupdate_args) +{ + // return immediately if no healty leds + if (!_overall_health) { + return; + } + + // get semaphore + _state_desired_semaphore = true; + + // check for all instances + if (paramupdate_args->instance == OREOLED_INSTANCE_ALL) { + // store desired pattern for all LEDs + for (uint8_t i = 0; i < OREOLED_NUM_LEDS; i++) { + if (_state_desired[i].mode != OREOLED_MODE_PATTERN_PARAM) { + _state_desired[i].mode = OREOLED_MODE_PATTERN_PARAM; + memcpy(&_desired_param_update[i], paramupdate_args, sizeof(_desired_param_update[0])); + _desired_param_update[i].instance = i; + } + } + _send_required = true; + } else if (paramupdate_args->instance < OREOLED_NUM_LEDS) { + // store desired pattern for one LED + if (_state_desired[paramupdate_args->instance].mode != OREOLED_MODE_PATTERN_PARAM) { + _state_desired[paramupdate_args->instance].mode = OREOLED_MODE_PATTERN_PARAM; + memcpy(&_desired_param_update[paramupdate_args->instance], paramupdate_args, sizeof(_desired_param_update[0])); + } + _send_required = true; + } + + // release semaphore + _state_desired_semaphore = false; +} + // set_rgb - set color as a combination of red, green and blue values for one or all LEDs void OreoLED_PX4::set_rgb(uint8_t instance, uint8_t red, uint8_t green, uint8_t blue) { @@ -334,7 +407,10 @@ void OreoLED_PX4::update_timer(void) if (!(_state_desired[i] == _state_sent[i])) { switch (_state_desired[i].mode) { case OREOLED_MODE_PATTERN: - // not yet supported + ioctl(_oreoled_fd, OREOLED_SET_PATTERN, (unsigned long)&_desired_pattern[i]); + break; + case OREOLED_MODE_PATTERN_PARAM: + ioctl(_oreoled_fd, OREOLED_UPDATE_PARAM, (unsigned long)&_desired_param_update[i]); break; case OREOLED_MODE_MACRO: { @@ -349,10 +425,13 @@ void OreoLED_PX4::update_timer(void) } break; case OREOLED_MODE_SYNC: - { ioctl(_oreoled_fd, OREOLED_FORCE_SYNC, 0); - } break; + default: + break; + } + if (_mavlink_override) { + _state_desired[i].mode = OREOLED_MODE_OVERRIDE; } // save state change _state_sent[i] = _state_desired[i]; @@ -371,29 +450,83 @@ void OreoLED_PX4::handle_led_control(mavlink_message_t *msg) return; } - // decode mavlink message - mavlink_led_control_t packet; - mavlink_msg_led_control_decode(msg, &packet); + _mavlink_override = true; - // exit immediately if instance is invalid - if (packet.instance >= OREOLED_NUM_LEDS && packet.instance != OREOLED_INSTANCE_ALL) { - return; - } + switch (msg->msgid) { + case MAVLINK_MSG_ID_LED_CONTROL_PATTERN: { + // decode mavlink message + mavlink_led_control_pattern_t packet; + mavlink_msg_led_control_pattern_decode(msg, &packet); - // if pattern is OFF, we clear pattern override so normal lighting should resume - if (packet.pattern == LED_CONTROL_PATTERN_OFF) { - _pattern_override = 0; - return; - } + // exit immediately if instance is invalid + if (packet.instance >= OREOLED_NUM_LEDS && packet.instance != OREOLED_INSTANCE_ALL) { + return; + } - // custom patterns not implemented - if (packet.pattern == LED_CONTROL_PATTERN_CUSTOM) { - return; - } + // handle the special "stop" pattern which returns LED control to AP_Notify + if (packet.pattern == LED_CONTROL_PATTERN_STOP) { + _mavlink_override = false; + return; + } + + // build the set pattern struct from the mavlink packet + oreoled_patternset_t setpattern; + setpattern.instance = packet.instance; + setpattern.pattern = (oreoled_pattern)packet.pattern; + setpattern.bias_red = packet.bias_red; + setpattern.bias_green = packet.bias_green; + setpattern.bias_blue = packet.bias_blue; + setpattern.amplitude_red = packet.amplitude_red; + setpattern.amplitude_green = packet.amplitude_green; + setpattern.amplitude_blue = packet.amplitude_blue; + setpattern.period = packet.period; + setpattern.repeat = packet.repeat; + setpattern.phase_offset = packet.phase_offset; + + set_pattern(&setpattern); + _mavlink_override = true; + } + break; + + case MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM: { + // decode mavlink message + mavlink_led_control_pattern_param_t packet; + mavlink_msg_led_control_pattern_param_decode(msg, &packet); + + // exit immediately if instance is invalid + if (packet.instance >= OREOLED_NUM_LEDS && packet.instance != OREOLED_INSTANCE_ALL) { + return; + } - // other patterns sent as macro - set_macro(packet.instance, (oreoled_macro)packet.pattern); - _pattern_override = packet.pattern; + // build the param update struct from the mavlink packet + oreoled_paramupdate_t paramupdate; + paramupdate.instance = packet.instance; + paramupdate.param = (oreoled_param)packet.param_type; + paramupdate.value = packet.param_value; + + set_pattern_param(¶mupdate); + _mavlink_override = true; + } + break; + + case MAVLINK_MSG_ID_LED_CONTROL_MACRO: { + // decode mavlink message + mavlink_led_control_macro_t packet; + mavlink_msg_led_control_macro_decode(msg, &packet); + + // exit immediately if instance is invalid + if (packet.instance >= OREOLED_NUM_LEDS && packet.instance != OREOLED_INSTANCE_ALL) { + return; + } + + set_macro(packet.instance, (oreoled_macro)packet.macro); + _mavlink_override = true; + } + break; + + default: + break; + } } #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_Notify/OreoLED_PX4.h b/libraries/AP_Notify/OreoLED_PX4.h index ff923a1cc9..d14ad94a5c 100644 --- a/libraries/AP_Notify/OreoLED_PX4.h +++ b/libraries/AP_Notify/OreoLED_PX4.h @@ -43,13 +43,19 @@ class OreoLED_PX4 : public NotifyDevice // healthy - return true if at least one LED is responding bool healthy() const { return _overall_health; } - // handle a LED_CONTROL message, by default device ignore message + // handle a LED_CONTROL messages void handle_led_control(mavlink_message_t *msg); private: // update_timer - called by scheduler and updates PX4 driver with commands void update_timer(void); + // set_pattern - set a pattern with all parameters + void set_pattern(oreoled_patternset_t *pattern_args); + + // set_pattern_param - set an individual pattern parameter + void set_pattern_param(oreoled_paramupdate_t *paramupdate_args); + // set_rgb - set color as a combination of red, green and blue values for one or all LEDs void set_rgb(uint8_t instance, uint8_t red, uint8_t green, uint8_t blue); @@ -59,9 +65,11 @@ class OreoLED_PX4 : public NotifyDevice // send_sync - force a syncronisation of the LEDs void send_sync(void); - // oreo led modes (pattern, macro or rgb) + // oreo led modes enum oreoled_mode { + OREOLED_MODE_OVERRIDE, OREOLED_MODE_PATTERN, + OREOLED_MODE_PATTERN_PARAM, OREOLED_MODE_MACRO, OREOLED_MODE_RGB, OREOLED_MODE_SYNC @@ -78,7 +86,8 @@ class OreoLED_PX4 : public NotifyDevice // operator== inline bool operator==(const oreo_state &os) { - return ((os.mode==mode) && (os.pattern==pattern) && (os.macro==macro) && (os.red==red) && (os.green==green) && (os.blue==blue)); + return ((os.mode==mode) && (os.pattern==pattern) && (os.macro==macro) && + (os.red==red) && (os.green==green) && (os.blue==blue)); } }; @@ -89,7 +98,9 @@ class OreoLED_PX4 : public NotifyDevice volatile bool _state_desired_semaphore; // true when we are updating the state desired values to ensure they are not sent prematurely oreo_state _state_desired[OREOLED_NUM_LEDS]; // desired state oreo_state _state_sent[OREOLED_NUM_LEDS]; // last state sent to led - uint8_t _pattern_override; // holds last processed pattern override, 0 if we are not overriding a pattern + oreoled_patternset_t _desired_pattern[OREOLED_NUM_LEDS]; + oreoled_paramupdate_t _desired_param_update[OREOLED_NUM_LEDS]; + bool _mavlink_override; // flag indicating if the LED is being overridden by mavlink }; #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index 9892c42c2c..2b1b486885 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -16,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 0, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 0, 0, 0, 0, 0, 0, 36, 60, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 40, 2, 206, 7, 29, 0, 0, 0, 0, 27, 44, 22, 0, 0, 0, 0, 0, 0, 42, 14, 2, 3, 2, 1, 33, 1, 6, 2, 4, 2, 3, 2, 8, 3, 3, 6, 7, 2, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 0, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 0, 0, 0, 0, 0, 0, 36, 60, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 40, 2, 206, 7, 15, 6, 4, 0, 0, 27, 44, 22, 0, 0, 0, 0, 0, 0, 42, 14, 2, 3, 2, 1, 33, 1, 6, 2, 4, 2, 3, 2, 8, 3, 3, 6, 7, 2, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 0, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 0, 0, 0, 0, 0, 0, 154, 178, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 229, 85, 159, 186, 72, 0, 0, 0, 0, 92, 36, 71, 0, 0, 0, 0, 0, 0, 134, 205, 94, 128, 54, 63, 112, 201, 221, 226, 238, 103, 235, 14, 69, 101, 50, 202, 17, 162, 0, 0, 0, 0, 0, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 0, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 0, 0, 0, 0, 0, 0, 154, 178, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 229, 85, 159, 186, 87, 101, 39, 0, 0, 92, 36, 71, 0, 0, 0, 0, 0, 0, 134, 205, 94, 128, 54, 63, 112, 201, 221, 226, 238, 103, 235, 14, 69, 101, 50, 202, 17, 162, 0, 0, 0, 0, 0, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"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_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, {"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_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"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_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, MAVLINK_MESSAGE_INFO_BATTERY2, MAVLINK_MESSAGE_INFO_AHRS3, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST, MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK, MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS, MAVLINK_MESSAGE_INFO_LED_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_MAG_CAL_PROGRESS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_GIMBAL_REPORT, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL, MAVLINK_MESSAGE_INFO_GIMBAL_RESET, MAVLINK_MESSAGE_INFO_GIMBAL_AXIS_CALIBRATION_PROGRESS, MAVLINK_MESSAGE_INFO_GIMBAL_SET_HOME_OFFSETS, MAVLINK_MESSAGE_INFO_GIMBAL_HOME_OFFSET_CALIBRATION_RESULT, MAVLINK_MESSAGE_INFO_GIMBAL_SET_FACTORY_PARAMETERS, MAVLINK_MESSAGE_INFO_GIMBAL_FACTORY_PARAMETERS_LOADED, MAVLINK_MESSAGE_INFO_GIMBAL_ERASE_FIRMWARE_AND_CONFIG, MAVLINK_MESSAGE_INFO_GIMBAL_PERFORM_FACTORY_TESTS, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT_FACTORY_TESTS_PROGRESS, MAVLINK_MESSAGE_INFO_GIMBAL_REQUEST_AXIS_CALIBRATION_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT_AXIS_CALIBRATION_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_REQUEST_AXIS_CALIBRATION, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT, MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT, MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE, MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_GPS_ACCURACY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"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_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, {"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_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"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_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, MAVLINK_MESSAGE_INFO_BATTERY2, MAVLINK_MESSAGE_INFO_AHRS3, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST, MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK, MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS, MAVLINK_MESSAGE_INFO_LED_CONTROL_PATTERN, MAVLINK_MESSAGE_INFO_LED_CONTROL_PATTERN_PARAM, MAVLINK_MESSAGE_INFO_LED_CONTROL_MACRO, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_GIMBAL_REPORT, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL, MAVLINK_MESSAGE_INFO_GIMBAL_RESET, MAVLINK_MESSAGE_INFO_GIMBAL_AXIS_CALIBRATION_PROGRESS, MAVLINK_MESSAGE_INFO_GIMBAL_SET_HOME_OFFSETS, MAVLINK_MESSAGE_INFO_GIMBAL_HOME_OFFSET_CALIBRATION_RESULT, MAVLINK_MESSAGE_INFO_GIMBAL_SET_FACTORY_PARAMETERS, MAVLINK_MESSAGE_INFO_GIMBAL_FACTORY_PARAMETERS_LOADED, MAVLINK_MESSAGE_INFO_GIMBAL_ERASE_FIRMWARE_AND_CONFIG, MAVLINK_MESSAGE_INFO_GIMBAL_PERFORM_FACTORY_TESTS, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT_FACTORY_TESTS_PROGRESS, MAVLINK_MESSAGE_INFO_GIMBAL_REQUEST_AXIS_CALIBRATION_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT_AXIS_CALIBRATION_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_REQUEST_AXIS_CALIBRATION, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT, MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT, MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE, MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_GPS_ACCURACY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -565,15 +565,69 @@ typedef enum GOPRO_BURST_RATE #endif /** @brief */ -#ifndef HAVE_ENUM_LED_CONTROL_PATTERN -#define HAVE_ENUM_LED_CONTROL_PATTERN -typedef enum LED_CONTROL_PATTERN +#ifndef HAVE_ENUM_LED_POSITIONS +#define HAVE_ENUM_LED_POSITIONS +typedef enum LED_POSITIONS { - LED_CONTROL_PATTERN_OFF=0, /* LED patterns off (return control to regular vehicle control) | */ - LED_CONTROL_PATTERN_FIRMWAREUPDATE=1, /* LEDs show pattern during firmware update | */ - LED_CONTROL_PATTERN_CUSTOM=255, /* Custom Pattern using custom bytes fields | */ - LED_CONTROL_PATTERN_ENUM_END=256, /* | */ -} LED_CONTROL_PATTERN; + LED_POSITION_BACK_LEFT=0, /* | */ + LED_POSITION_BACK_RIGHT=1, /* | */ + LED_POSITION_FRONT_RIGHT=2, /* | */ + LED_POSITION_FRONT_LEFT=3, /* | */ + LED_POSITION_ALL=255, /* | */ + LED_POSITIONS_ENUM_END=256, /* | */ +} LED_POSITIONS; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_LED_CONTROL_PATTERNS +#define HAVE_ENUM_LED_CONTROL_PATTERNS +typedef enum LED_CONTROL_PATTERNS +{ + LED_CONTROL_PATTERN_OFF=0, /* | */ + LED_CONTROL_PATTERN_BREATHE=1, /* | */ + LED_CONTROL_PATTERN_SOLID=2, /* | */ + LED_CONTROL_PATTERN_SIREN=3, /* | */ + LED_CONTROL_PATTERN_STROBE=4, /* | */ + LED_CONTROL_PATTERN_AVIATION_STROBE=5, /* | */ + LED_CONTROL_PATTERN_FADEIN=6, /* | */ + LED_CONTROL_PATTERN_FADEOUT=7, /* | */ + LED_CONTROL_PATTERN_STOP=255, /* LED patterns off (return control to regular vehicle control) | */ + LED_CONTROL_PATTERNS_ENUM_END=256, /* | */ +} LED_CONTROL_PATTERNS; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_LED_CONTROL_PARAMS +#define HAVE_ENUM_LED_CONTROL_PARAMS +typedef enum LED_CONTROL_PARAMS +{ + LED_CONTROL_PARAM_BIAS_RED=0, /* Bias of the red LED brightness | */ + LED_CONTROL_PARAM_BIAS_GREEN=1, /* Bias of the green LED brightness | */ + LED_CONTROL_PARAM_BIAS_BLUE=2, /* Bias of the blue LED brightness | */ + LED_CONTROL_PARAM_AMPLITUDE_RED=3, /* Amplitude of the red LED brightness | */ + LED_CONTROL_PARAM_AMPLITUDE_GREEN=4, /* Amplitude of the green LED brightness | */ + LED_CONTROL_PARAM_AMPLITUDE_BLUE=5, /* Amplitude of the blue LED brightness | */ + LED_CONTROL_PARAM_PERIOD=6, /* Pattern period (milliseconds) | */ + LED_CONTROL_PARAM_REPEAT=7, /* Numer of pattern cycles to run | */ + LED_CONTROL_PARAM_PHASEOFFSET=8, /* Pattern phase-offset (degrees) | */ + LED_CONTROL_PARAMS_ENUM_END=9, /* | */ +} LED_CONTROL_PARAMS; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_LED_CONTROL_MACROS +#define HAVE_ENUM_LED_CONTROL_MACROS +typedef enum LED_CONTROL_MACROS +{ + LED_CONTROL_MACRO_FWUPDATE=1, /* | */ + LED_CONTROL_MACRO_BREATHE=2, /* | */ + LED_CONTROL_MACRO_FADE_OUT=3, /* | */ + LED_CONTROL_MACRO_AMBER=4, /* | */ + LED_CONTROL_MACRO_WHITE=5, /* | */ + LED_CONTROL_MACRO_AUTOMOBILE=6, /* | */ + LED_CONTROL_MACRO_AVIATION=7, /* | */ + LED_CONTROL_MACROS_ENUM_END=8, /* | */ +} LED_CONTROL_MACROS; #endif /** @brief Flags in EKF_STATUS message */ @@ -681,7 +735,9 @@ typedef enum MAV_REMOTE_LOG_DATA_BLOCK_STATUSES #include "./mavlink_msg_autopilot_version_request.h" #include "./mavlink_msg_remote_log_data_block.h" #include "./mavlink_msg_remote_log_block_status.h" -#include "./mavlink_msg_led_control.h" +#include "./mavlink_msg_led_control_pattern.h" +#include "./mavlink_msg_led_control_pattern_param.h" +#include "./mavlink_msg_led_control_macro.h" #include "./mavlink_msg_mag_cal_progress.h" #include "./mavlink_msg_mag_cal_report.h" #include "./mavlink_msg_ekf_status_report.h" diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control.h deleted file mode 100644 index 42f7c1f2c7..0000000000 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control.h +++ /dev/null @@ -1,321 +0,0 @@ -// MESSAGE LED_CONTROL PACKING - -#define MAVLINK_MSG_ID_LED_CONTROL 186 - -typedef struct __mavlink_led_control_t -{ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t instance; /*< Instance (LED instance to control or 255 for all LEDs)*/ - uint8_t pattern; /*< Pattern (see LED_PATTERN_ENUM)*/ - uint8_t custom_len; /*< Custom Byte Length*/ - uint8_t custom_bytes[24]; /*< Custom Bytes*/ -} mavlink_led_control_t; - -#define MAVLINK_MSG_ID_LED_CONTROL_LEN 29 -#define MAVLINK_MSG_ID_186_LEN 29 - -#define MAVLINK_MSG_ID_LED_CONTROL_CRC 72 -#define MAVLINK_MSG_ID_186_CRC 72 - -#define MAVLINK_MSG_LED_CONTROL_FIELD_CUSTOM_BYTES_LEN 24 - -#define MAVLINK_MESSAGE_INFO_LED_CONTROL { \ - "LED_CONTROL", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_t, target_component) }, \ - { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_t, instance) }, \ - { "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_t, pattern) }, \ - { "custom_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_t, custom_len) }, \ - { "custom_bytes", NULL, MAVLINK_TYPE_UINT8_T, 24, 5, offsetof(mavlink_led_control_t, custom_bytes) }, \ - } \ -} - - -/** - * @brief Pack a led_control 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 target_system System ID - * @param target_component Component ID - * @param instance Instance (LED instance to control or 255 for all LEDs) - * @param pattern Pattern (see LED_PATTERN_ENUM) - * @param custom_len Custom Byte Length - * @param custom_bytes Custom Bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_led_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, instance); - _mav_put_uint8_t(buf, 3, pattern); - _mav_put_uint8_t(buf, 4, custom_len); - _mav_put_uint8_t_array(buf, 5, custom_bytes, 24); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#else - mavlink_led_control_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.instance = instance; - packet.pattern = pattern; - packet.custom_len = custom_len; - mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LED_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a led_control 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 target_system System ID - * @param target_component Component ID - * @param instance Instance (LED instance to control or 255 for all LEDs) - * @param pattern Pattern (see LED_PATTERN_ENUM) - * @param custom_len Custom Byte Length - * @param custom_bytes Custom Bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_led_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t instance,uint8_t pattern,uint8_t custom_len,const uint8_t *custom_bytes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, instance); - _mav_put_uint8_t(buf, 3, pattern); - _mav_put_uint8_t(buf, 4, custom_len); - _mav_put_uint8_t_array(buf, 5, custom_bytes, 24); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#else - mavlink_led_control_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.instance = instance; - packet.pattern = pattern; - packet.custom_len = custom_len; - mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LED_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a led_control 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 led_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_led_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_t* led_control) -{ - return mavlink_msg_led_control_pack(system_id, component_id, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes); -} - -/** - * @brief Encode a led_control 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 led_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_led_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_t* led_control) -{ - return mavlink_msg_led_control_pack_chan(system_id, component_id, chan, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes); -} - -/** - * @brief Send a led_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param instance Instance (LED instance to control or 255 for all LEDs) - * @param pattern Pattern (see LED_PATTERN_ENUM) - * @param custom_len Custom Byte Length - * @param custom_bytes Custom Bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_led_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, instance); - _mav_put_uint8_t(buf, 3, pattern); - _mav_put_uint8_t(buf, 4, custom_len); - _mav_put_uint8_t_array(buf, 5, custom_bytes, 24); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -#else - mavlink_led_control_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.instance = instance; - packet.pattern = pattern; - packet.custom_len = custom_len; - mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LED_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient 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_led_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, instance); - _mav_put_uint8_t(buf, 3, pattern); - _mav_put_uint8_t(buf, 4, custom_len); - _mav_put_uint8_t_array(buf, 5, custom_bytes, 24); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -#else - mavlink_led_control_t *packet = (mavlink_led_control_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->instance = instance; - packet->pattern = pattern; - packet->custom_len = custom_len; - mav_array_memcpy(packet->custom_bytes, custom_bytes, sizeof(uint8_t)*24); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LED_CONTROL UNPACKING - - -/** - * @brief Get field target_system from led_control message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_led_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from led_control message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_led_control_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field instance from led_control message - * - * @return Instance (LED instance to control or 255 for all LEDs) - */ -static inline uint8_t mavlink_msg_led_control_get_instance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field pattern from led_control message - * - * @return Pattern (see LED_PATTERN_ENUM) - */ -static inline uint8_t mavlink_msg_led_control_get_pattern(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field custom_len from led_control message - * - * @return Custom Byte Length - */ -static inline uint8_t mavlink_msg_led_control_get_custom_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field custom_bytes from led_control message - * - * @return Custom Bytes - */ -static inline uint16_t mavlink_msg_led_control_get_custom_bytes(const mavlink_message_t* msg, uint8_t *custom_bytes) -{ - return _MAV_RETURN_uint8_t_array(msg, custom_bytes, 24, 5); -} - -/** - * @brief Decode a led_control message into a struct - * - * @param msg The message to decode - * @param led_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_led_control_decode(const mavlink_message_t* msg, mavlink_led_control_t* led_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - led_control->target_system = mavlink_msg_led_control_get_target_system(msg); - led_control->target_component = mavlink_msg_led_control_get_target_component(msg); - led_control->instance = mavlink_msg_led_control_get_instance(msg); - led_control->pattern = mavlink_msg_led_control_get_pattern(msg); - led_control->custom_len = mavlink_msg_led_control_get_custom_len(msg); - mavlink_msg_led_control_get_custom_bytes(msg, led_control->custom_bytes); -#else - memcpy(led_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LED_CONTROL_LEN); -#endif -} diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_macro.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_macro.h new file mode 100644 index 0000000000..457b83325f --- /dev/null +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_macro.h @@ -0,0 +1,281 @@ +// MESSAGE LED_CONTROL_MACRO PACKING + +#define MAVLINK_MSG_ID_LED_CONTROL_MACRO 188 + +typedef struct __mavlink_led_control_macro_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t instance; /*< Instance (see LED_POSITIONS)*/ + uint8_t macro; /*< Pattern (see LED_CONTROL_MACROS)*/ +} mavlink_led_control_macro_t; + +#define MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN 4 +#define MAVLINK_MSG_ID_188_LEN 4 + +#define MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC 39 +#define MAVLINK_MSG_ID_188_CRC 39 + + + +#define MAVLINK_MESSAGE_INFO_LED_CONTROL_MACRO { \ + "LED_CONTROL_MACRO", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_macro_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_macro_t, target_component) }, \ + { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_macro_t, instance) }, \ + { "macro", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_macro_t, macro) }, \ + } \ +} + + +/** + * @brief Pack a led_control_macro 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param macro Pattern (see LED_CONTROL_MACROS) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_macro_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t macro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, instance); + _mav_put_uint8_t(buf, 3, macro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#else + mavlink_led_control_macro_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.macro = macro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_MACRO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +} + +/** + * @brief Pack a led_control_macro 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param macro Pattern (see LED_CONTROL_MACROS) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_macro_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t instance,uint8_t macro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, instance); + _mav_put_uint8_t(buf, 3, macro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#else + mavlink_led_control_macro_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.macro = macro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_MACRO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +} + +/** + * @brief Encode a led_control_macro 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 led_control_macro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_macro_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_macro_t* led_control_macro) +{ + return mavlink_msg_led_control_macro_pack(system_id, component_id, msg, led_control_macro->target_system, led_control_macro->target_component, led_control_macro->instance, led_control_macro->macro); +} + +/** + * @brief Encode a led_control_macro 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 led_control_macro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_macro_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_macro_t* led_control_macro) +{ + return mavlink_msg_led_control_macro_pack_chan(system_id, component_id, chan, msg, led_control_macro->target_system, led_control_macro->target_component, led_control_macro->instance, led_control_macro->macro); +} + +/** + * @brief Send a led_control_macro message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param macro Pattern (see LED_CONTROL_MACROS) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_led_control_macro_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t macro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, instance); + _mav_put_uint8_t(buf, 3, macro); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +#else + mavlink_led_control_macro_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.macro = macro; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient 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_led_control_macro_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t macro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, instance); + _mav_put_uint8_t(buf, 3, macro); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, buf, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +#else + mavlink_led_control_macro_t *packet = (mavlink_led_control_macro_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + packet->instance = instance; + packet->macro = macro; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN, MAVLINK_MSG_ID_LED_CONTROL_MACRO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_MACRO, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LED_CONTROL_MACRO UNPACKING + + +/** + * @brief Get field target_system from led_control_macro message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_led_control_macro_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from led_control_macro message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_led_control_macro_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field instance from led_control_macro message + * + * @return Instance (see LED_POSITIONS) + */ +static inline uint8_t mavlink_msg_led_control_macro_get_instance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field macro from led_control_macro message + * + * @return Pattern (see LED_CONTROL_MACROS) + */ +static inline uint8_t mavlink_msg_led_control_macro_get_macro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a led_control_macro message into a struct + * + * @param msg The message to decode + * @param led_control_macro C-struct to decode the message contents into + */ +static inline void mavlink_msg_led_control_macro_decode(const mavlink_message_t* msg, mavlink_led_control_macro_t* led_control_macro) +{ +#if MAVLINK_NEED_BYTE_SWAP + led_control_macro->target_system = mavlink_msg_led_control_macro_get_target_system(msg); + led_control_macro->target_component = mavlink_msg_led_control_macro_get_target_component(msg); + led_control_macro->instance = mavlink_msg_led_control_macro_get_instance(msg); + led_control_macro->macro = mavlink_msg_led_control_macro_get_macro(msg); +#else + memcpy(led_control_macro, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LED_CONTROL_MACRO_LEN); +#endif +} diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern.h new file mode 100644 index 0000000000..da7edaf634 --- /dev/null +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern.h @@ -0,0 +1,497 @@ +// MESSAGE LED_CONTROL_PATTERN PACKING + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN 186 + +typedef struct __mavlink_led_control_pattern_t +{ + uint16_t period; /*< Pattern period (milliseconds)*/ + uint16_t phase_offset; /*< Pattern phase-offset (degrees)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t instance; /*< Instance (see LED_POSITIONS)*/ + uint8_t pattern; /*< Pattern (see LED_CONTROL_PATTERNS)*/ + uint8_t bias_red; /*< Bias of the red LED brightness*/ + uint8_t bias_green; /*< Bias of the green LED brightness*/ + uint8_t bias_blue; /*< Bias of the blue LED brightness*/ + uint8_t amplitude_red; /*< Amplitude of the red LED brightness*/ + uint8_t amplitude_green; /*< Amplitude of the green LED brightness*/ + uint8_t amplitude_blue; /*< Amplitude of the blue LED brightness*/ + int8_t repeat; /*< Numer of pattern cycles to run*/ +} mavlink_led_control_pattern_t; + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN 15 +#define MAVLINK_MSG_ID_186_LEN 15 + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC 87 +#define MAVLINK_MSG_ID_186_CRC 87 + + + +#define MAVLINK_MESSAGE_INFO_LED_CONTROL_PATTERN { \ + "LED_CONTROL_PATTERN", \ + 13, \ + { { "period", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_led_control_pattern_t, period) }, \ + { "phase_offset", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_led_control_pattern_t, phase_offset) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_pattern_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_led_control_pattern_t, target_component) }, \ + { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_led_control_pattern_t, instance) }, \ + { "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_led_control_pattern_t, pattern) }, \ + { "bias_red", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_led_control_pattern_t, bias_red) }, \ + { "bias_green", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_led_control_pattern_t, bias_green) }, \ + { "bias_blue", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_led_control_pattern_t, bias_blue) }, \ + { "amplitude_red", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_led_control_pattern_t, amplitude_red) }, \ + { "amplitude_green", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_led_control_pattern_t, amplitude_green) }, \ + { "amplitude_blue", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_led_control_pattern_t, amplitude_blue) }, \ + { "repeat", NULL, MAVLINK_TYPE_INT8_T, 0, 14, offsetof(mavlink_led_control_pattern_t, repeat) }, \ + } \ +} + + +/** + * @brief Pack a led_control_pattern 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param pattern Pattern (see LED_CONTROL_PATTERNS) + * @param bias_red Bias of the red LED brightness + * @param bias_green Bias of the green LED brightness + * @param bias_blue Bias of the blue LED brightness + * @param amplitude_red Amplitude of the red LED brightness + * @param amplitude_green Amplitude of the green LED brightness + * @param amplitude_blue Amplitude of the blue LED brightness + * @param period Pattern period (milliseconds) + * @param repeat Numer of pattern cycles to run + * @param phase_offset Pattern phase-offset (degrees) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_pattern_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t bias_red, uint8_t bias_green, uint8_t bias_blue, uint8_t amplitude_red, uint8_t amplitude_green, uint8_t amplitude_blue, uint16_t period, int8_t repeat, uint16_t phase_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN]; + _mav_put_uint16_t(buf, 0, period); + _mav_put_uint16_t(buf, 2, phase_offset); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, instance); + _mav_put_uint8_t(buf, 7, pattern); + _mav_put_uint8_t(buf, 8, bias_red); + _mav_put_uint8_t(buf, 9, bias_green); + _mav_put_uint8_t(buf, 10, bias_blue); + _mav_put_uint8_t(buf, 11, amplitude_red); + _mav_put_uint8_t(buf, 12, amplitude_green); + _mav_put_uint8_t(buf, 13, amplitude_blue); + _mav_put_int8_t(buf, 14, repeat); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#else + mavlink_led_control_pattern_t packet; + packet.period = period; + packet.phase_offset = phase_offset; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.pattern = pattern; + packet.bias_red = bias_red; + packet.bias_green = bias_green; + packet.bias_blue = bias_blue; + packet.amplitude_red = amplitude_red; + packet.amplitude_green = amplitude_green; + packet.amplitude_blue = amplitude_blue; + packet.repeat = repeat; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_PATTERN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +} + +/** + * @brief Pack a led_control_pattern 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param pattern Pattern (see LED_CONTROL_PATTERNS) + * @param bias_red Bias of the red LED brightness + * @param bias_green Bias of the green LED brightness + * @param bias_blue Bias of the blue LED brightness + * @param amplitude_red Amplitude of the red LED brightness + * @param amplitude_green Amplitude of the green LED brightness + * @param amplitude_blue Amplitude of the blue LED brightness + * @param period Pattern period (milliseconds) + * @param repeat Numer of pattern cycles to run + * @param phase_offset Pattern phase-offset (degrees) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_pattern_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t instance,uint8_t pattern,uint8_t bias_red,uint8_t bias_green,uint8_t bias_blue,uint8_t amplitude_red,uint8_t amplitude_green,uint8_t amplitude_blue,uint16_t period,int8_t repeat,uint16_t phase_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN]; + _mav_put_uint16_t(buf, 0, period); + _mav_put_uint16_t(buf, 2, phase_offset); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, instance); + _mav_put_uint8_t(buf, 7, pattern); + _mav_put_uint8_t(buf, 8, bias_red); + _mav_put_uint8_t(buf, 9, bias_green); + _mav_put_uint8_t(buf, 10, bias_blue); + _mav_put_uint8_t(buf, 11, amplitude_red); + _mav_put_uint8_t(buf, 12, amplitude_green); + _mav_put_uint8_t(buf, 13, amplitude_blue); + _mav_put_int8_t(buf, 14, repeat); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#else + mavlink_led_control_pattern_t packet; + packet.period = period; + packet.phase_offset = phase_offset; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.pattern = pattern; + packet.bias_red = bias_red; + packet.bias_green = bias_green; + packet.bias_blue = bias_blue; + packet.amplitude_red = amplitude_red; + packet.amplitude_green = amplitude_green; + packet.amplitude_blue = amplitude_blue; + packet.repeat = repeat; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_PATTERN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +} + +/** + * @brief Encode a led_control_pattern 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 led_control_pattern C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_pattern_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_pattern_t* led_control_pattern) +{ + return mavlink_msg_led_control_pattern_pack(system_id, component_id, msg, led_control_pattern->target_system, led_control_pattern->target_component, led_control_pattern->instance, led_control_pattern->pattern, led_control_pattern->bias_red, led_control_pattern->bias_green, led_control_pattern->bias_blue, led_control_pattern->amplitude_red, led_control_pattern->amplitude_green, led_control_pattern->amplitude_blue, led_control_pattern->period, led_control_pattern->repeat, led_control_pattern->phase_offset); +} + +/** + * @brief Encode a led_control_pattern 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 led_control_pattern C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_pattern_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_pattern_t* led_control_pattern) +{ + return mavlink_msg_led_control_pattern_pack_chan(system_id, component_id, chan, msg, led_control_pattern->target_system, led_control_pattern->target_component, led_control_pattern->instance, led_control_pattern->pattern, led_control_pattern->bias_red, led_control_pattern->bias_green, led_control_pattern->bias_blue, led_control_pattern->amplitude_red, led_control_pattern->amplitude_green, led_control_pattern->amplitude_blue, led_control_pattern->period, led_control_pattern->repeat, led_control_pattern->phase_offset); +} + +/** + * @brief Send a led_control_pattern message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param pattern Pattern (see LED_CONTROL_PATTERNS) + * @param bias_red Bias of the red LED brightness + * @param bias_green Bias of the green LED brightness + * @param bias_blue Bias of the blue LED brightness + * @param amplitude_red Amplitude of the red LED brightness + * @param amplitude_green Amplitude of the green LED brightness + * @param amplitude_blue Amplitude of the blue LED brightness + * @param period Pattern period (milliseconds) + * @param repeat Numer of pattern cycles to run + * @param phase_offset Pattern phase-offset (degrees) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_led_control_pattern_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t bias_red, uint8_t bias_green, uint8_t bias_blue, uint8_t amplitude_red, uint8_t amplitude_green, uint8_t amplitude_blue, uint16_t period, int8_t repeat, uint16_t phase_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN]; + _mav_put_uint16_t(buf, 0, period); + _mav_put_uint16_t(buf, 2, phase_offset); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, instance); + _mav_put_uint8_t(buf, 7, pattern); + _mav_put_uint8_t(buf, 8, bias_red); + _mav_put_uint8_t(buf, 9, bias_green); + _mav_put_uint8_t(buf, 10, bias_blue); + _mav_put_uint8_t(buf, 11, amplitude_red); + _mav_put_uint8_t(buf, 12, amplitude_green); + _mav_put_uint8_t(buf, 13, amplitude_blue); + _mav_put_int8_t(buf, 14, repeat); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +#else + mavlink_led_control_pattern_t packet; + packet.period = period; + packet.phase_offset = phase_offset; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.pattern = pattern; + packet.bias_red = bias_red; + packet.bias_green = bias_green; + packet.bias_blue = bias_blue; + packet.amplitude_red = amplitude_red; + packet.amplitude_green = amplitude_green; + packet.amplitude_blue = amplitude_blue; + packet.repeat = repeat; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient 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_led_control_pattern_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t bias_red, uint8_t bias_green, uint8_t bias_blue, uint8_t amplitude_red, uint8_t amplitude_green, uint8_t amplitude_blue, uint16_t period, int8_t repeat, uint16_t phase_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, period); + _mav_put_uint16_t(buf, 2, phase_offset); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, instance); + _mav_put_uint8_t(buf, 7, pattern); + _mav_put_uint8_t(buf, 8, bias_red); + _mav_put_uint8_t(buf, 9, bias_green); + _mav_put_uint8_t(buf, 10, bias_blue); + _mav_put_uint8_t(buf, 11, amplitude_red); + _mav_put_uint8_t(buf, 12, amplitude_green); + _mav_put_uint8_t(buf, 13, amplitude_blue); + _mav_put_int8_t(buf, 14, repeat); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +#else + mavlink_led_control_pattern_t *packet = (mavlink_led_control_pattern_t *)msgbuf; + packet->period = period; + packet->phase_offset = phase_offset; + packet->target_system = target_system; + packet->target_component = target_component; + packet->instance = instance; + packet->pattern = pattern; + packet->bias_red = bias_red; + packet->bias_green = bias_green; + packet->bias_blue = bias_blue; + packet->amplitude_red = amplitude_red; + packet->amplitude_green = amplitude_green; + packet->amplitude_blue = amplitude_blue; + packet->repeat = repeat; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LED_CONTROL_PATTERN UNPACKING + + +/** + * @brief Get field target_system from led_control_pattern message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from led_control_pattern message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field instance from led_control_pattern message + * + * @return Instance (see LED_POSITIONS) + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_instance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field pattern from led_control_pattern message + * + * @return Pattern (see LED_CONTROL_PATTERNS) + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_pattern(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field bias_red from led_control_pattern message + * + * @return Bias of the red LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_bias_red(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field bias_green from led_control_pattern message + * + * @return Bias of the green LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_bias_green(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field bias_blue from led_control_pattern message + * + * @return Bias of the blue LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_bias_blue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field amplitude_red from led_control_pattern message + * + * @return Amplitude of the red LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_amplitude_red(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field amplitude_green from led_control_pattern message + * + * @return Amplitude of the green LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_amplitude_green(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field amplitude_blue from led_control_pattern message + * + * @return Amplitude of the blue LED brightness + */ +static inline uint8_t mavlink_msg_led_control_pattern_get_amplitude_blue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Get field period from led_control_pattern message + * + * @return Pattern period (milliseconds) + */ +static inline uint16_t mavlink_msg_led_control_pattern_get_period(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field repeat from led_control_pattern message + * + * @return Numer of pattern cycles to run + */ +static inline int8_t mavlink_msg_led_control_pattern_get_repeat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 14); +} + +/** + * @brief Get field phase_offset from led_control_pattern message + * + * @return Pattern phase-offset (degrees) + */ +static inline uint16_t mavlink_msg_led_control_pattern_get_phase_offset(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a led_control_pattern message into a struct + * + * @param msg The message to decode + * @param led_control_pattern C-struct to decode the message contents into + */ +static inline void mavlink_msg_led_control_pattern_decode(const mavlink_message_t* msg, mavlink_led_control_pattern_t* led_control_pattern) +{ +#if MAVLINK_NEED_BYTE_SWAP + led_control_pattern->period = mavlink_msg_led_control_pattern_get_period(msg); + led_control_pattern->phase_offset = mavlink_msg_led_control_pattern_get_phase_offset(msg); + led_control_pattern->target_system = mavlink_msg_led_control_pattern_get_target_system(msg); + led_control_pattern->target_component = mavlink_msg_led_control_pattern_get_target_component(msg); + led_control_pattern->instance = mavlink_msg_led_control_pattern_get_instance(msg); + led_control_pattern->pattern = mavlink_msg_led_control_pattern_get_pattern(msg); + led_control_pattern->bias_red = mavlink_msg_led_control_pattern_get_bias_red(msg); + led_control_pattern->bias_green = mavlink_msg_led_control_pattern_get_bias_green(msg); + led_control_pattern->bias_blue = mavlink_msg_led_control_pattern_get_bias_blue(msg); + led_control_pattern->amplitude_red = mavlink_msg_led_control_pattern_get_amplitude_red(msg); + led_control_pattern->amplitude_green = mavlink_msg_led_control_pattern_get_amplitude_green(msg); + led_control_pattern->amplitude_blue = mavlink_msg_led_control_pattern_get_amplitude_blue(msg); + led_control_pattern->repeat = mavlink_msg_led_control_pattern_get_repeat(msg); +#else + memcpy(led_control_pattern, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LED_CONTROL_PATTERN_LEN); +#endif +} diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern_param.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern_param.h new file mode 100644 index 0000000000..be7fc965fd --- /dev/null +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_led_control_pattern_param.h @@ -0,0 +1,305 @@ +// MESSAGE LED_CONTROL_PATTERN_PARAM PACKING + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM 187 + +typedef struct __mavlink_led_control_pattern_param_t +{ + uint16_t param_value; /*< Parameter value*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t instance; /*< Instance (see LED_POSITIONS)*/ + uint8_t param_type; /*< Parameter type (see LED_CONTROL_PARAMS)*/ +} mavlink_led_control_pattern_param_t; + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN 6 +#define MAVLINK_MSG_ID_187_LEN 6 + +#define MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC 101 +#define MAVLINK_MSG_ID_187_CRC 101 + + + +#define MAVLINK_MESSAGE_INFO_LED_CONTROL_PATTERN_PARAM { \ + "LED_CONTROL_PATTERN_PARAM", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_led_control_pattern_param_t, param_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_pattern_param_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_pattern_param_t, target_component) }, \ + { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_pattern_param_t, instance) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_led_control_pattern_param_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a led_control_pattern_param 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param param_type Parameter type (see LED_CONTROL_PARAMS) + * @param param_value Parameter value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_pattern_param_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t param_type, uint16_t param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN]; + _mav_put_uint16_t(buf, 0, param_value); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, instance); + _mav_put_uint8_t(buf, 5, param_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#else + mavlink_led_control_pattern_param_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.param_type = param_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +} + +/** + * @brief Pack a led_control_pattern_param 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 target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param param_type Parameter type (see LED_CONTROL_PARAMS) + * @param param_value Parameter value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_led_control_pattern_param_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t instance,uint8_t param_type,uint16_t param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN]; + _mav_put_uint16_t(buf, 0, param_value); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, instance); + _mav_put_uint8_t(buf, 5, param_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#else + mavlink_led_control_pattern_param_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.param_type = param_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +} + +/** + * @brief Encode a led_control_pattern_param 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 led_control_pattern_param C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_pattern_param_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_pattern_param_t* led_control_pattern_param) +{ + return mavlink_msg_led_control_pattern_param_pack(system_id, component_id, msg, led_control_pattern_param->target_system, led_control_pattern_param->target_component, led_control_pattern_param->instance, led_control_pattern_param->param_type, led_control_pattern_param->param_value); +} + +/** + * @brief Encode a led_control_pattern_param 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 led_control_pattern_param C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_led_control_pattern_param_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_pattern_param_t* led_control_pattern_param) +{ + return mavlink_msg_led_control_pattern_param_pack_chan(system_id, component_id, chan, msg, led_control_pattern_param->target_system, led_control_pattern_param->target_component, led_control_pattern_param->instance, led_control_pattern_param->param_type, led_control_pattern_param->param_value); +} + +/** + * @brief Send a led_control_pattern_param message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param instance Instance (see LED_POSITIONS) + * @param param_type Parameter type (see LED_CONTROL_PARAMS) + * @param param_value Parameter value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_led_control_pattern_param_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t param_type, uint16_t param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN]; + _mav_put_uint16_t(buf, 0, param_value); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, instance); + _mav_put_uint8_t(buf, 5, param_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +#else + mavlink_led_control_pattern_param_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.instance = instance; + packet.param_type = param_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient 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_led_control_pattern_param_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t param_type, uint16_t param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, param_value); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, instance); + _mav_put_uint8_t(buf, 5, param_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, buf, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +#else + mavlink_led_control_pattern_param_t *packet = (mavlink_led_control_pattern_param_t *)msgbuf; + packet->param_value = param_value; + packet->target_system = target_system; + packet->target_component = target_component; + packet->instance = instance; + packet->param_type = param_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LED_CONTROL_PATTERN_PARAM UNPACKING + + +/** + * @brief Get field target_system from led_control_pattern_param message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_led_control_pattern_param_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from led_control_pattern_param message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_led_control_pattern_param_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field instance from led_control_pattern_param message + * + * @return Instance (see LED_POSITIONS) + */ +static inline uint8_t mavlink_msg_led_control_pattern_param_get_instance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field param_type from led_control_pattern_param message + * + * @return Parameter type (see LED_CONTROL_PARAMS) + */ +static inline uint8_t mavlink_msg_led_control_pattern_param_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_value from led_control_pattern_param message + * + * @return Parameter value + */ +static inline uint16_t mavlink_msg_led_control_pattern_param_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a led_control_pattern_param message into a struct + * + * @param msg The message to decode + * @param led_control_pattern_param C-struct to decode the message contents into + */ +static inline void mavlink_msg_led_control_pattern_param_decode(const mavlink_message_t* msg, mavlink_led_control_pattern_param_t* led_control_pattern_param) +{ +#if MAVLINK_NEED_BYTE_SWAP + led_control_pattern_param->param_value = mavlink_msg_led_control_pattern_param_get_param_value(msg); + led_control_pattern_param->target_system = mavlink_msg_led_control_pattern_param_get_target_system(msg); + led_control_pattern_param->target_component = mavlink_msg_led_control_pattern_param_get_target_component(msg); + led_control_pattern_param->instance = mavlink_msg_led_control_pattern_param_get_instance(msg); + led_control_pattern_param->param_type = mavlink_msg_led_control_pattern_param_get_param_type(msg); +#else + memcpy(led_control_pattern_param, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LED_CONTROL_PATTERN_PARAM_LEN); +#endif +} diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 785313fee1..e59ac623a4 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -1704,38 +1704,45 @@ static void mavlink_test_remote_log_block_status(uint8_t system_id, uint8_t comp MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } -static void mavlink_test_led_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +static void mavlink_test_led_control_pattern(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) { mavlink_message_t msg; uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; - mavlink_led_control_t packet_in = { - 5,72,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107 } + mavlink_led_control_pattern_t packet_in = { + 17235,17339,17,84,151,218,29,96,163,230,41,108,175 }; - mavlink_led_control_t packet1, packet2; + mavlink_led_control_pattern_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); + packet1.period = packet_in.period; + packet1.phase_offset = packet_in.phase_offset; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; packet1.instance = packet_in.instance; packet1.pattern = packet_in.pattern; - packet1.custom_len = packet_in.custom_len; + packet1.bias_red = packet_in.bias_red; + packet1.bias_green = packet_in.bias_green; + packet1.bias_blue = packet_in.bias_blue; + packet1.amplitude_red = packet_in.amplitude_red; + packet1.amplitude_green = packet_in.amplitude_green; + packet1.amplitude_blue = packet_in.amplitude_blue; + packet1.repeat = packet_in.repeat; - mav_array_memcpy(packet1.custom_bytes, packet_in.custom_bytes, sizeof(uint8_t)*24); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_led_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_led_control_decode(&msg, &packet2); + mavlink_msg_led_control_pattern_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_led_control_pattern_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_led_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.custom_len , packet1.custom_bytes ); - mavlink_msg_led_control_decode(&msg, &packet2); + mavlink_msg_led_control_pattern_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.bias_red , packet1.bias_green , packet1.bias_blue , packet1.amplitude_red , packet1.amplitude_green , packet1.amplitude_blue , packet1.period , packet1.repeat , packet1.phase_offset ); + mavlink_msg_led_control_pattern_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_led_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.custom_len , packet1.custom_bytes ); - mavlink_msg_led_control_decode(&msg, &packet2); + mavlink_msg_led_control_pattern_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.bias_red , packet1.bias_green , packet1.bias_blue , packet1.amplitude_red , packet1.amplitude_green , packet1.amplitude_blue , packet1.period , packet1.repeat , packet1.phase_offset ); + mavlink_msg_led_control_pattern_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); @@ -1743,12 +1750,105 @@ static void mavlink_test_led_control(uint8_t system_id, uint8_t component_id, ma for (i=0; i - - - LED patterns off (return control to regular vehicle control) - LEDs show pattern during firmware update - Custom Pattern using custom bytes fields + + + + + + + + + + + + + + + + + + + + + LED patterns off (return control to regular vehicle control) + + + + + + + Bias of the red LED brightness + + + Bias of the green LED brightness + + + Bias of the blue LED brightness + + + Amplitude of the red LED brightness + + + Amplitude of the green LED brightness + + + Amplitude of the blue LED brightness + + + Pattern period (milliseconds) + + + Numer of pattern cycles to run + + + Pattern phase-offset (degrees) + + + + + + + + + + + + @@ -1152,14 +1211,38 @@ log data block status - - Control vehicle LEDs + + Control vehicle LED brightness pattern + System ID + Component ID + Instance (see LED_POSITIONS) + Pattern (see LED_CONTROL_PATTERNS) + Bias of the red LED brightness + Bias of the green LED brightness + Bias of the blue LED brightness + Amplitude of the red LED brightness + Amplitude of the green LED brightness + Amplitude of the blue LED brightness + Pattern period (milliseconds) + Numer of pattern cycles to run + Pattern phase-offset (degrees) + + + + Control vehicle LED pattern parameters + System ID + Component ID + Instance (see LED_POSITIONS) + Parameter type (see LED_CONTROL_PARAMS) + Parameter value + + + + Control vehicle LED predefined macros System ID Component ID - Instance (LED instance to control or 255 for all LEDs) - Pattern (see LED_PATTERN_ENUM) - Custom Byte Length - Custom Bytes + Instance (see LED_POSITIONS) + Pattern (see LED_CONTROL_MACROS) diff --git a/mk/PX4/ROMFS/firmware/oreoled.bin b/mk/PX4/ROMFS/firmware/oreoled.bin index a8b058b2e8..b6e52d8bb1 100644 Binary files a/mk/PX4/ROMFS/firmware/oreoled.bin and b/mk/PX4/ROMFS/firmware/oreoled.bin differ